Note: This tutorial refers to software in the electric distribution.. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Planning Description Configuration Wizard
Description: This tutorial explains the use of the planning description configuration wizard, which automatically generates a stack containing configuration and launch files used in arm planning.Keywords: planning, wizard, ros, arm, navigation, electric
Tutorial Level: INTERMEDIATE
Next Tutorial: Understanding the Autogenerated Arm Navigation Application Planning Components Visualizer
Introduction
One of the primary goals of the 1.0 release of arm navigation in E-Turtle is to make it easier to use the software on new manipulators. To that end we have developed a tool that creates an arm navigation application given a URDF description file. Towards this end we have developed a wizard application - the Planning Description Configuration Wizard - that will guide you through the creation of your arm navigation application.
At the end of this tutorial you will have done the following for your robot:
- Set up the planning groups - primarily kinematic chains for manipulators - for your robot.
- Generated the setup for testing for self-collisions of robot links
- Generated launch files for numerical inverse kinematics solvers for your kinematic chain
- Generated configuration for randomized joint space planners and trajectory filters for your planning groups
- Generated launch files for an application that will allow to view the different components of the arm navigation system and an application that should actually execute collision-free trajectories when attached to your mechanism controllers.
Prerequisites
The primary prerequisite for this tutorial is that you have a URDF file for your robot. In order to create this file you should follow one of the URDF tutorials. Once you have a URDF file for your robot, make sure that it is fully expanded from the .xacro format to the .xml format. If the resulting file does not have a warning like the following you probably haven't done the conversion correctly:
<!-- ==================================================================== --> <!-- | This document was autogenerated by xacro from pr2.urdf.xacro | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- =================================================================-->
Your URDF file should exist in a ros package in the $ROS_PACKAGE_PATH of your system, and all of your resources (including meshes and materials) should be available in this package. The wizard will use the collision models (added under the <collision> tag in the URDF) if they are available. Otherwise it will use the <visual> tag geometry.
You also must have installed the package 'ros-electric-arm-navigation' and its prerequisites.
You can run this tutorial for the PR2 by using test files contained in the arm navigation stack in the package planning_models directory test_urdf. We will be using this as an example throughout this tutorial.
Launching The Wizard
Attention: As this will load Rviz with a new configuration, be sure to have saved your old config. You might even rescue it from ~/.rviz/ if the 'bad' Rviz is still running.
To launch the wizard, open up a terminal and enter the following:
roslaunch planning_environment planning_description_configuration_wizard.launch urdf_package:=<Your urdf package name> urdf_path:=<relative path to the urdf file in your urdf package>
This will bring up an Rviz window with the proper configuration, and a window containing the wizard itself. In Rviz, you should see your robot's visual URDF model and a planar grid. The wizard is designed to run alongside Rviz, and interacting with the wizard will display markers in Rviz.
To run the wizard with the PR2 use the following command:
roslaunch planning_environment planning_description_configuration_wizard.launch urdf_package:=planning_models urdf_path:=test_urdf/robot.xml
Using The Wizard
The wizard is a graphical program which should guide you through the automatic generation of a set of configuration and launch files for your robot. The first step of the wizard is to choose a configuration mode, and a sampling mode.
The Initial Configuration Screen
There are two decisions you must make on the initial screen of the wizard. For most users "Easy" mode and the "Normal" setting for sampling density should be used.
Configuration Modes
The wizard has two modes: an "Easy" mode, and an "Advanced" mode. In "Easy" mode, the wizard will automatically generate configuration files without much intervention on your part, while the "Advanced" mode allows you to manually configure a number of different parts of the configuration process. If it's your first time using the wizard use the easy mode.
Sampling Modes
To generate configuration files for your robot, the wizard will automatically sample a large number of joint states, and check the robot for self collisions in these states. With more samples, the wizard can generate a more accurate picture of your robot's kinematic properties. The wizard provides five sampling densities, from "Very Dense" to "Very Sparse." To get the most accurate results you can use a denser sampling, but the program can take a very long time to run (on the order of hours). Sparser sampling methods will go very quickly, from minutes down to seconds.
Planning Groups (Easy and Advanced Mode)
In either mode the most important part of the configuration is creating your planning groups. Planning groups are groupings of parts of your robot that you are interested in using in arm navigation applications. For instance, if you have a single arm on your robot with a manipulator on the end that arm will need its own planning group.
Once you've selected a configuration mode and a sampling mode, you can move on to selecting planning groups by pressing "Next". The wizard provides two methods of creating planning groups: Kinematic Chains and Joint Collections. To access these methods press either the "Add Kinematic Chain Group" button or the "Add Joint Collection Group" button. You must have at least one valid group to proceed through the wizard - if you don't have a valid group the "Done with groups" button at the bottom will be greyed out. Note that most robots will only have kinematic chain groups - one for each manipulator. Arm navigation may have trouble generating plans for arbitrary joint collections.
Kinematic Chains
A kinematic chain for a robot is a series of joints and links in your robot tree that follow a direct path of ancestry. For our purposes a kinematic chain is configured by a selecting a base link and a tip link. The kinematic chain is determined by starting at the tip link and traversing up the kinematic tree until the base link is reached - the traversed joints and links make up the planning group. For a manipulator the tip link of a kinematic chain is typically the end effector link (excluding grippers or fingers) of the robot, while the base link is typically a link fixed to the base of the robot. If the base link cannot be reached by traversing up the kinematic tree from the tip link then the kinematic chain is not valid.
In the planning group selection window, you will see a tree representing all of the links in your robot and their connections to one another. By clicking the arrows next to names you can expand further levels of the tree. You can also just type link names directly into the text boxes if you already know what they should be. When you select a link in the tree the corresponding link should be highlighted with blue lines in Rviz. Select the base link, and tip link from this tree structure, name your planning group, and press the "Add Group" button. The wizard will validate your new planning group to ensure that it is a valid kinematic chain. If the group is valid it will appear as markers in Rviz. Verify that all the links of your chain are colored green and that the end effector is colored in magenta. Warning you may need to set an alpha value lower than 1.0 in your robot model to see the link colors. At this point you can return to the group menu, stay on this page, or advance to the next stage of the configuration process. If you get informed that there's an error be sure that you are setting your base and tip links such that they represent a valid kinematic chain and try to add the group again.
For the PR2 we configured the right arm as shown:
And Rviz shows the following (with a lower alpha in the robot model):
Joint Collections
A joint collection is an arbitrary group of joints that form a planning group for the robot. Inverse kinematics is not necessarily defined for a group of joints, and we will not configure IK for these groups, but the planning can still potentially plan in joint space for them.
At the joint collections page, you can select an arbitrary group of joints to be in your planning group. Your group must be named and consist of at least one link - once you have done with you can add the group using the "Add Group" button. The links that are part of the joint collection will be shown in Rviz in green, and all links lower on the kinematic tree will be shown in magenta.
After adding a joint collection group you will have the option to remain on this page, return to the group page, or proceed with the configuration.
Advanced Mode options
These options are only available in advanced mode - most users won't need to use them.
A Note on Determining Self-collision Operations
One of the primary things this program does is to attempt to determine which pairs of links in your robot's body should have collision checking enabled or disabled during self-collision checking. Self-collision checking is very important - generating plans that cause the robot to collide with itself can result in damage to the robot. Our randomized planners depend on having reliable binary self-collision checking during the search for a motion plan - they must be able to test whether a configuration results in harmful collision between different links of the robot. One of the complicating factors is that some parts of the robot's body can naturally and safely be in collision with each other - any two links that meet at a joint will likely geometrically intersect without causing issues.
Our system functions by first assuming that all collisions are harmful. We then determine the pairs of links that need not be checked for collision. There are two classes of link pairs for which we would like to disable collisions. The first and most important are link pairs that are always or frequently in collision by design, but can collide safely. Links that are adjacent or near each other in the robot and will always or frequently be in collision belong to this group. We need to disable these collision pairs to get accurate binary collision checking - if we detect self-collision in all or virtually all states our planners will not be able to function. Our secondary goal is to make self-collision checking as fast as possible - the bulk of the computation cost of determining a plan is determining whether or not states are in collision, so we would like to reduce the time required for doing this check. Thus we would also like to distinguish pairs of links that can never be in collision with each other - where collision is physically impossible. This is especially important for situations where link pairs are physically near each other but can't contact. In these cases if we fail to disable collision checking for this pair then every time we test for self-collision we will need to do a costly collision test for those pairs; this takes time and is unnecessary for safety.
The method we use to try to determine which link pairs belong to these two classes is to sample randomly in the full joint space of your robot - picking random values in the legal joint limits for each joint - and then get the full list of colliding link pairs for each resulting state. We then track the incidence of collision between links and attempt to classify different link pairs: whether links are adjacent, are always or frequently in collision, whether they are in collision in the default state, and whether they are never in collision. In the advanced mode we allow you to change the behavior of the sampling and provide options to change the default behavior.
Degree of Freedom Selection
If you are running the wizard in advanced mode, then after selecting planning groups, the wizard will prompt you to select degrees of freedom to sample during the collision checking process. Enabled joints will be run through their limits during collision checking, while disabled joints will remain in their default states. By default all joints are enabled. Even advanced users will not generally need to alter these values.
Reducing the number of joints sampled during the self-collision classification process will help focus on the parts of the joint space that affect collisions most. For instance, your robot may have high-degree of freedom hands that you aren't planning to directly motion plan for. By disabling those joints for sampling you will leave them in the default state, and the search space will be narrowed to include only those joints which are important to sample. Additionally, if you have a number of joints in the base of your robot that will not affect self-collisions then these joints can be safely disabled. On the PR2 all of the caster joints fall under this categorization.
Adjacent Links
The next screen you will encounter in advanced mode will show you all the adjacent links in your robot's kinematic tree. Links that are separated by a single joint are said to be adjacent. By default self-collision checking between these link pairs is disabled, but in advanced mode these collisions can be selectively enabled. If you have two adjacent links that should be tested for self-collision enable that collision check here. If you elect to disable adjacent pairs that link pair will not be considered in future tests.
Other Self Collision Categories
The next several screens walk you through the process of categorization of different kinds of collision pairs. First we determine links that are always in collision - these links are found to be in collision in every sampled pose. These collisions are disabled - arm navigation will not be able to function with them enabled.
We next check for collisions when the robot is in the default joint state. The default state. The default state for a single-DOF joint is specified as 0.0 if that is a valid value for the joint - otherwise, the default value is the midpoint between the lower and upper joint limits. You can optionally enable or disable these collisions.
We next look for pairs that are in collision a high percentage of the time - in 50% or more of the samples. Having such high incidence of self-collision is going to make it more time consuming to plan for your robot. These link pairs are disabled by default.
The final classification is the most time consuming - in this test we attempt to distinguish between link pairs that cannot possibly be in collision and those that can be in collision even if the incidence is very rare. The more dense the sampling the more accurate the differentiation between these two classes. The output for this stage will be lists of pairs that collide and those that don't, with collision incidence rates for those pairs that do collide. Clicking on a colliding pair will show the pose and the site of the pairwise collision in Rviz. You can customize which pairs will and will not be checked for collisions - by default any link pairs that collide in any samples will be enabled by default, and pairs that never collide will have collision checking disabled.
Wizard file output
In either Easy or Advanced mode you will finally be prompted for a location to put your new application package - note that a full ROS package will be created, and it's most convenient to select a location within a stack that's already in your ROS package path so that you can get access to your application easily. The package name will be "<your_robot_name>_arm_navigation." Note that the program will remove any directory of the same name in your chosen parent directory. Note that you must make sure that your preferred parent location or the individual package location are included in the $ROS_PACKAGE_PATH environment variable.
For more information on the contents of your new application, as well as things in the application you may want to configure, see the tutorial on Understanding the Autogenerated Arm Navigation Application.
To start visually experimenting with the components that arm navigation makes available for your robot see the tutorial on the Planning Components Visualizer